Skip to content


ardupilot  None  ros2  dds  micro ros  xrce  lua  sitl  scripts  plugin  gazebo  garden  SITL  debug  rangefinder  pymavlink  mavros  distance sensor  system_time  timesync  ardurover  script  cheat sheet  mavlink  wireshark  mavproxy  mission planner  cmake  gtest  ctest  101  cpp  c++  format  fmt  smart pointers  multithreading  spdlog  cyclonedds  eprosima  fastdds  aptly  apt  repository  repo  local  mirror  encryption  pgp  docker  arm  container  state  networking  network  nvidia  python  app  devcontainer  gui  tutorial  tips  volume  mount  compose  multi-stage  stage  docker compose  microsoft  dotnet  .net  c#  vscode  git  bundle  backup  submodules  github  hooks  pre-commit  marpit  presentation  marp  markdown  mermaid  mkdocs  qml  qt  qtcreator  video  ffmpeg  gstreamer  cheat-sheet  sdp  opencv  appsrc  appsink  acceleration  va-api  intel  v4l2loopback  pipe  compositor  alpha  shmsink  shmsrc  intersink  intersrc  tee  queue  udp  stream  gst  binding  gi  kml  geo  gis  spatial  gdal  ogr  raster  vector  qgc  qgroundcontrol  snippets  cheat Sheet  asyncio  event  future  thread  task  can  canbus  click  cli  cupy  numpy  gpu  dataclass  slots  dev container  fastapi  rest  uvicorn  deb  debian  package  setup  stdeb  project  jupyter  widgets  interactive  plot  matplotlib  ipywidgets  3d  subplot  open3d  point cloud  template  black  isort  templates  cookiecutter  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  from a-z  fixture  scope  logging  pytest.ini  mock  parameterize  enum  flag  iterator  generator  yaml  yml  logging config  tuple  namedtuple  typing  annotation  generic  literal  protocol  self  typed dict  typevar  pyzmq  zmq  msgpack  slam  cartographer  slam_toolbox  action  namespace  remap  control2  demo  diff-drive  ignition  ros2_control  effort  velocity  gdb  qos  tag  plugins  msg  node  zero-copy  shm  rmw  discovery  zenoh  bridge  zenoh-plugin-ros2dds  algorithm  calibration  diff  pid  dev  colcon  colcon_cd  clean  custom  bloom  settings  behavior  py_trees  bt  behavior_trees  blackboard  visualization  debugging  diagnostic  DiagnosticTask  diagnostics  tutorials  math  apm  rat_runtime_monitor  bag  rosbag  rosbags  tools  ros  smach  state machine  web  rosbridge  vue  profile  gazebo-classic  launch  spawn  model  cook  camera  sensors  gps  imu  ray  gazebo_ros_ray_sensor  lidar  ultrsonic  range  ultrasonic  gazebo classic  wrench  gazebo_ros_state  gz  sdf  world  vscode tips  gazebogz-sim-joint-position-controller-system  simulation  ros_gz_bridge  ign  xacro  diff_drive  odom  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  tmuxp  nav  nav2  turtlebot  perception  test  rclpy  goal abort  cancel goal  action client  action server  custom messages  executor  MultiThreadedExecutor  SingleThreadedExecutor  lifecycle  parameter  param  dynamic-reconfigure  get  global server  persist_parameter  service  client  setup.py  package.xml  parameters  msgs  executers  pub  sub  rqt  rviz  rviz2  pose  marker  tf2  local_setup  rosdep  package manager  project settings  vcstool  urdf  robot_state_publisher  urdf_to_graphiz  joint  link  rust  deep learning  ai  beginner  regression  reinforcement learning  q learning  gym  gymnasium  deepsort  onnx  inference  build  source  wheel  cuda  vision  siam-mask  tracking  segmentation  yolo  ultralytics  yolov8  jetson  tensorrt  rest api  js  javascript  async  cross-compiler  esp32  nano  i2c  adafruit  arduino  sensor  mb1202  uart  serial  tfmini  gpio  embedded  rpi  raspberry pi  arducam  teensy  microros  udev  rule  usb  micro python  pymakr  config  material  workshope  texture  joints  loop device  rootfs  zah  linux  rm  ubuntu  sudo  sudoers  nopasswd  visudo  shell  key  gpg  sign  commands  update-alternative  dpkg  ip  ss  netstat  snap  deploy  ssh  systemd  socat  tc  mtu  select  robotics  path planning  trajectory  speed  pcl  kalman_filter  kalman  filter  control  code  extensions  remote  json  schema  yocto  poky  qemu  projects  courses to follow  matrix  graphics  rotation  2d  course  drone  quad  uav  geometric control  se3  so3  joint_states  JointState  Header  vrx  buoyancy 

Part8 - QoS

ROS2 QoS allows users to fine-tune the transmission behavior according to their own applications


Topics in ROS2 have three dimensions:

  • Name: string
  • Type: msg type like std_msgs/String
  • QoS: Define extra promises about the pub/sub behavior

QoS#

  • QoS Policy: QoS “type” or “setting”
  • QoS Profile: A complete group of all policies
  • QoS Offer:
  • QoS Request:
  • Compatibility:
check topic qos settings
ros2 topic info --verbose </topic name>

Policy#

Policy Description
History Keep last: only store up to N samples, configurable via the queue depth option.
Keep all: store all samples, subject to the configured resource limits of the underlying middleware.
Depth Depth of history queue when specifying Keep last
Reliability Best effort: attempt to deliver samples, but may lose them if the network is not robust.
Reliable: guarantee that samples are delivered, may retry multiple times.
Durability Transient local: the publisher becomes responsible for persisting samples for “late-joining” subscribers.
Volatile: no attempt is made to persist samples.
Deadline Duration: the expected maximum amount of time between subsequent messages being published to a topic
Lifespan how long the sent message can live
Liveliness Liveliness sets the Lease Duration, and the publisher is considered offline after a certain time
Automatic
Manual by topic

Profile#

A QoS profile defines a set of policies that are expected to go well together for a particular use case.
for example:

  • service_default
  • sensor_data
  • parameters
  • system_default

more info check ROS2 document

Sensor data#

For sensor data, in most cases it’s more important to receive readings in a timely fashion, rather than ensuring that all of them arrive. That is, developers want the latest samples as soon as they are captured, at the expense of maybe losing some. For that reason the sensor data profile uses best effort reliability and a smaller queue size.

profile define rmw_qos_profile_t

sensor_data
static const rmw_qos_profile_t rmw_qos_profile_sensor_data =
{
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
5,
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false
};

fields list

  • history
  • depth
  • reliability
  • durability
  • deadline
  • lifespan
  • liveliness
  • liveliness_lease_duration
  • avoid_ros_namespace_conventions

doc

Demos#

sub code pub cli#

  • Subscriber Node defined with sensor data QoS
  • Pub cli to publish message with compatibility QoS
subscriber
import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from std_msgs.msg import String

class MinimalSubQoS(Node):
    def __init__(self) -> None:
        super().__init__("minimal_sub_qos")

        self.__sub = self.create_subscription(
            String,
            "topic",
            self.__cb,
            qos_profile_sensor_data
        )
        self.__sub

    def __cb(self, msg:String):
        self.get_logger().info(msg.data)


def main(args=None):
    rclpy.init(args=args)
    sub_node = MinimalSubQoS()
    rclpy.spin(sub_node)
    sub_node.destroy_node()
    rclpy.shutdown()
pub cli
ros2 topic pub -1 --qos-profile sensor_data /topic std_msgs/msg/String "data: hello"

pub code sub cli#

publisher
import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from std_msgs.msg import String

class MinimalPubQos(Node):
    def __init__(self) -> None:
        super().__init__("minimal_pub_qos")

        self.__pub = self.create_publisher(
            String,
            "topic",
            qos_profile_sensor_data
        )
        self.__timer = self.create_timer(
            timer_period_sec=0.5,
            callback=self.__timer_cb)
        self.__counter = 0

    def __timer_cb(self):
        msg = String()
        msg.data = "Hello QoS {}".format(self.__counter)
        self.__pub.publish(msg)
        self.__counter += 1

def main(args=None):
    rclpy.init(args=args)
    pub_node = MinimalPubQos()
    rclpy.spin(pub_node)
    pub_node.destroy_node()
    rclpy.shutdown()
cli echo topic
# work
ros2 topic echo --qos-profile sensor_data /topic

# work
ros2 topic echo  /topic

# not work
ros2 topic echo --qos-profile services_default /topic

# work
ros2 topic echo --qos-reliability best_effort /topic

QoS compatibility#

In order for Publisher and Subscriber to establish a connection, the QoS set by the two must be compatible. DDS adopts the Request-Offer model. In short, the communication level provided by Publisher must be greater than or equal to that required by Subscriber. For detailed compatibility table, please refer to ROS2 official document


Reference#